Skip to content


ai  101  pytorch  classification  nvidia  cuda  install  tensorrt  yolo  ardupilot  None  ros2  dds  micro ros  xrce  sitl  plugin  SITL  debug  rangefinder  pymavlink  mavros  gazebo  distance sensor  system_time  timesync  cmake  gtest  ctest  cpp  c++  format  fmt  multithreading  spdlog  camera  coordinate system  orb  matching  opencv  build  transformation  computer vision  homography  optical flow  of  trackers  cv  cyclonedds  eprosima  fastdds  simulation  config  ignition  bridge  sdf  tips  ign-transport  sensors  lidar  aptly  apt  encryption  pgp  docker  git  bundle  github  hooks  pre-commit  lxd  container  lxc  x11  profile  vscode  marpit  presentation  marp  markdown  mermaid  video  ffmpeg  gstreamer  cheat-sheet  sdp  v4l2loopback  gi  snippets  cheat Sheet  python  asyncio  future  click  cli  numpy  project  template  black  isort  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  mock  iterator  generator  logging  tuple  namedtuple  typing  annotation  pyzmq  zmq  msgpack  action  namespace  remap  control2  ros2_control  gdb  qos  tag  plugins  msg  node  zero-copy  shm  tutorial  algorithm  calibration  diff  pid  dev  colcon  colcon_cd  rpi  arm  qemu  settings  behavior  plot  visualization  debugging  diagnostic  diagnostics  tutorials  gst  math  apm  rat_runtime_monitor  web  rosbridge  vue  binding  discovery  gazebo-classic  launch  spawn  cook  gps  imu  ray  gazebo_ros_ray_sensor  ultrsonic  range  ultrasonic  gazebo classic  wrench  effort  odom  ign  gz  xacro  ros_ign  diff_drive  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  nav  slam  test  rclpy  executor  MultiThreadedExecutor  SingleThreadedExecutor  param  dynamic-reconfigure  service  client  setup.py  package.xml  parameter  parameters  custom  msgs  executers  pub  sub  rqt  rviz  rviz2  pose  marker  tf2  deb  package  setup  local_setup  rosdep  package manager  project settings  vcstool  cross-compiler  nano  texture  tmuxp  rootfs  embedded  zah  linux  rm  ubuntu  ip  ss  network  netstat  snap  deploy  ssh  systemd  mkdocs  extensions  socat  networking  serial  udp  tc  mtu  select  px4  robotics  kalman_filter  kalman  filter  control  todo  vscode-ext  json  yaml  schema  yocto  poky  world  gazebo_ros2_control  position_controller  effort_controller  velocity_controller  urdf  gazebo_ros_force  gazebo_ros_joint_state_publisher  robot_state_publisher  joint_state_publisher  projects  vrx  buoyancy 

ROS2 rclpy executor#

By default, rclpy offers two different executors for the user to choose from:

  • SingleThreadedExecutor (default)
  • MultiThreadedExecutor

SingleThreadedExecutor: executes callbacks in a single thread, one at a time, and thus the previous callback must always finish before a new one can begin execution.

MultiThreadedExecutor: executing several callbacks simultaneously.

Callback groups#

ROS 2 allows organizing the callbacks of a node in groups.

  • MutuallyExclusiveCallbackGroup
  • ReentrantCallbackGroup

MutuallyExclusiveCallbackGroup: Callbacks of this group must not be executed in parallel.

ReentrantCallbackGroup: Callbacks of this group may be executed in parallel.

callback examples - subscription callback - timer callback - service callback (request on server) - action server and client callback - Future done callback

demo#

Node with timer that handle long time work, the demo assign timer callback to each type of group with MultiThreadedExecutor

ReentrantCallbackGroup#

ReentrantCallbackGroup
import rclpy
from rclpy.node import Node
from rclpy.executors import MultiThreadedExecutor
from rclpy.callback_groups import ReentrantCallbackGroup
import time
import threading

WORKER_THREAD = 10
WORKER_10HZ = 1/10
PAYLOAD_TIME = 1/2

class MyNode(Node):
    def __init__(self):
        node_name="executer_demo"
        super().__init__(node_name)
        g = ReentrantCallbackGroup()
        self.create_timer(WORKER_10HZ, self.__timer_handler, callback_group=g)
        self.get_logger().info("Hello ROS2")

    def __timer_handler(self):
        self.get_logger().info(f"work: {threading.current_thread().name}")
        time.sleep(PAYLOAD_TIME)

def main(args=None):
    rclpy.init(args=args)
    node = MyNode()
    try:
        exec = MultiThreadedExecutor(WORKER_THREAD)
        exec.add_node(node)
        exec.spin()
    except KeyboardInterrupt:
        print("User exit")
    finally:
        node.destroy_node()
        rclpy.try_shutdown()

if __name__ == '__main__':
    main()
[INFO] [1680619887.064644971] [keyboard]: work: ThreadPoolExecutor-0_2
[INFO] [1680619887.163538444] [keyboard]: work: ThreadPoolExecutor-0_3
[INFO] [1680619887.264196196] [keyboard]: work: ThreadPoolExecutor-0_4
[INFO] [1680619887.364816744] [keyboard]: work: ThreadPoolExecutor-0_5
[INFO] [1680619887.464378506] [keyboard]: work: ThreadPoolExecutor-0_0
[INFO] [1680619887.564040306] [keyboard]: work: ThreadPoolExecutor-0_6
[INFO] [1680619887.665020484] [keyboard]: work: ThreadPoolExecutor-0_1
[INFO] [1680619887.764469847] [keyboard]: work: ThreadPoolExecutor-0_2
[INFO] [1680619887.864734746] [keyboard]: work: ThreadPoolExecutor-0_3
[INFO] [1680619887.964096619] [keyboard]: work: ThreadPoolExecutor-0_4

The executer success to run payload in time interval 10hz

MutuallyExclusiveCallbackGroup#

MutuallyExclusiveCallbackGroup
import rclpy
from rclpy.node import Node
from rclpy.executors import MultiThreadedExecutor
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
import time
import threading

WORKER_THREAD = 10
WORKER_10HZ = 1/10
PAYLOAD_TIME = 1/2

class MyNode(Node):
    def __init__(self):
        node_name="executer_demo"
        super().__init__(node_name)
        g = MutuallyExclusiveCallbackGroup()
        self.create_timer(WORKER_10HZ, self.__timer_handler, callback_group=g)
        self.get_logger().info("Hello ROS2")

    def __timer_handler(self):
        self.get_logger().info(f"work: {threading.current_thread().name}")
        time.sleep(PAYLOAD_TIME)

def main(args=None):
    rclpy.init(args=args)
    node = MyNode()
    try:
        exec = MultiThreadedExecutor(WORKER_THREAD)
        exec.add_node(node)
        exec.spin()
    except KeyboardInterrupt:
        print("User exit")
    finally:
        node.destroy_node()
        rclpy.try_shutdown()

if __name__ == '__main__':
    main()
[INFO] [1680619992.063696171] [executer_demo]: work: ThreadPoolExecutor-0_0
[INFO] [1680619992.565431058] [executer_demo]: work: ThreadPoolExecutor-0_1
[INFO] [1680619993.068422713] [executer_demo]: work: ThreadPoolExecutor-0_0
[INFO] [1680619993.571697147] [executer_demo]: work: ThreadPoolExecutor-0_1
[INFO] [1680619994.073350571] [executer_demo]: work: ThreadPoolExecutor-0_0
[INFO] [1680619994.576600477] [executer_demo]: work: ThreadPoolExecutor-0_1

The timer success to run the payload only in serial one ofter anther#

Reference#